being.can package

All things CAN / CANopen.

Quick primer on CanOpen. CanOpen is a communication protocol that builds on top of CAN. There are two main ways of communication: SDO and PDO. The addresses for values are stored in the Object Dictionary with an index value and optionally with a sub-index. The index is commonly noted in hex.

There are many different standardized communication parameters device profiles. For motors of main interest are: - CiA 301 - CANopen application layer and communication profile - CiA 402 - CANopen device profile for drives and motion control

CiA 301 are some standard addresses. CiA 402 defines a device state machine, different operation modes, homing and communication procedure for triggering motion on the motors.

STORE_EDS: int = 0x1021

Some manufacturer use this for downloading the object dictionary directly from the device.

SUPPORTED_DEVICE_TYPES: Dict[bytes, str] = {b'\x92\x01\x02\x00': 'eds_files/maxon_EPOS4_50-5.eds', b'\x92\x01B\x00': 'eds_files/MCLM3002P-CO.eds'}

Device type bytes to local EDS file mapping.

sdo_client(network: canopen.network.Network, nodeId: int, od: Optional[canopen.objectdictionary.ObjectDictionary] = None) Iterator[canopen.sdo.client.SdoClient][source]

Temporary SDO client connection. Can be used for SDO communication connection without having an object dictionary / EDS at hand. Without object dictionary only integer based addresses are supported.

Parameters
  • network – Connected CANopen network.

  • nodeId – Node ID.

  • od (optional) – Object dictionary.

Yields

SdoClient instance.

Example

>>> with sdo_client(network, nodeId=8) as client:
...     deviceType = client.upload(0x1000, subindex=0)
load_object_dictionary(network: canopen.network.Network, nodeId: int) canopen.objectdictionary.ObjectDictionary[source]

Get object dictionary for node. Ping node, try to download EDS from it, see if we have a fallback. RuntimeError otherwise.

Parameters
  • network (Network / CanBackend) – Connected CAN network.

  • nodeId – Node ID to load object dictionary for.

Returns

Object dictionary for node.

Submodules

being.can.cia_301 module

CiA 301 object dictionary address definitions.

DEVICE_TYPE: int = 0x1000

Indication of the device type.

ERROR_REGISTER: int = 0x1001

Error register.

IDENTITY_OBJECT: int = 0x1018

Identity object.

VENDOR_ID: int = 1

Identity object vendor id subindex.

PRODUCT_CODE: int = 2

Identity object product code subindex.

REVISION_NUMBER: int = 3

Identity object revision number subindex.

SERIAL_NUMBER: int = 4

Identity object serial number subindex.

COB_ID_EMCY: int = 0x1014

CAN object identifier of the emergency object.

COB_ID_SYNC: int = 0x1005

CAN object identifier of the SYNC object.

MANUFACTURER_DEVICE_NAME: int = 0x1008

Device name.

MANUFACTURER_HARDWARE_VERSION: int = 0x1009

Hardware version.

MANUFACTURER_SOFTWARE_VERSION: int = 0x100a

Software version.

being.can.cia_402 module

CiA 402 object dictionary addresses, definitions, state machine and CiA402Node class.

CiA402Node is a trimmed down version of canopen.BaseNode402. We favor SDO communication during setup but synchronous acyclic PDO communication during operation. Also added support for being.can.cia_402.OperationMode.CYCLIC_SYNCHRONOUS_POSITION.

CONTROLWORD: int = 0x6040

Controlword.

STATUSWORD: int = 0x6041

Statusword.

MODES_OF_OPERATION: int = 0x6060

Selecting the active drive profile.

MODES_OF_OPERATION_DISPLAY: int = 0x6061

Get supported modes of operations for drive.

POSITION_DEMAND_VALUE: int = 0x6062

Target position in user units.

POSITION_ACTUAL_VALUE: int = 0x6064

Actual position in internal units.

POSITION_WINDOW: int = 0x6067

Target corridor around set-point value for target reached.

POSITION_WINDOW_TIME: int = 0x6068

Time needed in target corridor for target reached.

VELOCITY_DEMAND_VALUE: int = 0x606b

Target velocity in user units.

VELOCITY_ACTUAL_VALUE: int = 0x606c

Actual velocity in internal units.

TARGET_POSITION: int = 0x607a

Target position in internal units.

POSITION_RANGE_LIMIT: int = 0x607b

Min / max position range limit.

SOFTWARE_POSITION_LIMIT: int = 0x607d

Min / max software position range limit.

MIN_POSITION_LIMIT: int = 1

Subindex for lower position range limit.

MAX_POSITION_LIMIT: int = 2

Subindex for upper position range limit.

MAX_PROFILE_VELOCITY: int = 0x607f

Maximum velocity. Units vendor dependent.

PROFILE_VELOCITY: int = 0x6081

Maximum velocity. Units vendor dependent.

PROFILE_ACCELERATION: int = 0x6083

Maximum acceleration.

PROFILE_DECELERATION: int = 0x6084

Maximum deceleration.

QUICK_STOP_DECELERATION: int = 0x6085

Quick stop deceleration.

HOMING_METHOD: int = 0x6098

Homing method number.

HOMING_SPEEDS: int = 0x6099

Speed values of homing.

Homing speed for switch searching.

Homing speed for zero search.

HOMING_ACCELERATION: int = 0x609a

Acceleration during homing.

DIGITAL_INPUTS: int = 0x60fd

Read state of digital inputs (read-only).

TARGET_VELOCITY: int = 0x60ff

Target velocity.

SUPPORTED_DRIVE_MODES: int = 0x6502

Supported operating modes for drive.

class State(value)[source]

Bases: enum.Enum

CANopen CiA 402 states.

START = 1
NOT_READY_TO_SWITCH_ON = 2
SWITCH_ON_DISABLED = 3
READY_TO_SWITCH_ON = 4
SWITCHED_ON = 5
OPERATION_ENABLED = 6
QUICK_STOP_ACTIVE = 7
FAULT_REACTION_ACTIVE = 8
FAULT = 9
HALT = 10
class CW(value)[source]

Bases: enum.IntEnum

Controlword bits.

SWITCH_ON = 0b1
ENABLE_VOLTAGE = 0b10
QUICK_STOP = 0b100
ENABLE_OPERATION = 0b1000
NEW_SET_POINT = 0b10000
START_HOMING_OPERATION = 0b10000
ENABLE_IP_MODE = 0b10000
CHANGE_SET_IMMEDIATELY = 0b100000
ABS_REL = 0b1000000
FAULT_RESET = 0b10000000
HALT = 0b100000000
class Command(value)[source]

Bases: enum.IntEnum

CANopen CiA 402 controlword commands for state transitions.

SHUT_DOWN = 0b110
SWITCH_ON = 0b111
DISABLE_VOLTAGE = 0b0
QUICK_STOP = 0b10
DISABLE_OPERATION = 0b111
ENABLE_OPERATION = 0b1111
FAULT_RESET = 0b10000000
class SW(value)[source]

Bases: enum.IntEnum

Statusword bits.

READY_TO_SWITCH_ON = 0b1
SWITCHED_ON = 0b10
OPERATION_ENABLED = 0b100
FAULT = 0b1000
VOLTAGE_ENABLED = 0b10000
QUICK_STOP = 0b100000
SWITCH_ON_DISABLED = 0b1000000
WARNING = 0b10000000
REMOTE = 0b1000000000
TARGET_REACHED = 0b10000000000
INTERNAL_LIMIT_ACTIVE = 0b100000000000
ACKNOWLEDGE = 0b1000000000000
HOMING_ATTAINED = 0b1000000000000
HOMING_ERROR = 0b10000000000000
DEVIATION_ERROR = 0b10000000000000
class OperationMode(value)[source]

Bases: enum.IntEnum

Modes of Operation (0x6060 / 0x6061).

NO_MODE = 0
PROFILE_POSITION = 1
VELOCITY = 2
PROFILE_VELOCITY = 3
PROFILE_TORQUE = 4
HOMING = 6
INTERPOLATED_POSITION = 7
CYCLIC_SYNCHRONOUS_POSITION = 8
CYCLIC_SYNCHRONOUS_VELOCITY = 9
CYCLIC_SYNCHRONOUS_TORQUE = 10
OPEN_LOOP_SCALAR_MODE = -1
OPEN_LOOP_VECTOR_MODE = -2
TRANSITION_COMMANDS: Dict[Tuple[being.can.cia_402.State, being.can.cia_402.State], being.can.cia_402.Command]

Possible state transitions edges and the corresponding controlword command.

POSSIBLE_TRANSITIONS: Dict[being.can.cia_402.State, Set[being.can.cia_402.State]] = defaultdict(<class 'set'>, {<State.SWITCH_ON_DISABLED: 3>: {<State.READY_TO_SWITCH_ON: 4>}, <State.SWITCHED_ON: 5>: {<State.OPERATION_ENABLED: 6>, <State.READY_TO_SWITCH_ON: 4>, <State.SWITCH_ON_DISABLED: 3>}, <State.OPERATION_ENABLED: 6>: {<State.SWITCHED_ON: 5>, <State.QUICK_STOP_ACTIVE: 7>, <State.READY_TO_SWITCH_ON: 4>, <State.SWITCH_ON_DISABLED: 3>}, <State.READY_TO_SWITCH_ON: 4>: {<State.SWITCHED_ON: 5>, <State.SWITCH_ON_DISABLED: 3>}, <State.QUICK_STOP_ACTIVE: 7>: {<State.SWITCH_ON_DISABLED: 3>, <State.OPERATION_ENABLED: 6>}, <State.FAULT: 9>: {<State.SWITCH_ON_DISABLED: 3>}, <State.START: 1>: {<State.NOT_READY_TO_SWITCH_ON: 2>}, <State.NOT_READY_TO_SWITCH_ON: 2>: {<State.SWITCH_ON_DISABLED: 3>}, <State.FAULT_REACTION_ACTIVE: 8>: {<State.FAULT: 9>}, <State.HALT: 10>: set()})

Reachable states from a given start state.

VALID_OP_MODE_CHANGE_STATES: Set[being.can.cia_402.State] = {<State.READY_TO_SWITCH_ON: 4>, <State.SWITCH_ON_DISABLED: 3>, <State.SWITCHED_ON: 5>}

Not every state support switching of operation mode.

STATUSWORD_2_STATE: List[Tuple[int, int, being.can.cia_402.State]]

Statusword bit masks for state loopkup.

which_state(statusword: int) being.can.cia_402.State[source]

Extract state from statusword number.

Parameters

statusword – Statusword number.

Returns

Current state.

Raises

ValueError – If no valid state was found.

supported_operation_modes(supportedDriveModes: int) Iterator[being.can.cia_402.OperationMode][source]

Which operation modes are supported? Extract information from value of SUPPORTED_DRIVE_MODES (0x6502).

Parameters

supportedDriveModes – Received value from 0x6502.

Yields

Supported drive operation modes for the node.

POSITIVE: float = 1.0

Positive homing direction.

RISING: float = 1.0

Rising home switch edge.

NEGATIVE: float = -1.0

Negative direction.

FALLING: float = -1.0

Falling home switch edge.

UNAVAILABLE: float = 0.0

Unavailable indicator.

UNDEFINED: float = 0.0

Undefined indicator.

class HomingParam(endSwitch: float = 0.0, homeSwitch: float = 0.0, homeSwitchEdge: float = 0.0, indexPulse: bool = False, direction: float = 0.0, hardStop: bool = False)[source]

Bases: NamedTuple

Intermediate homing parameters representation to describe the different CiA 402 homing methods.

Create new instance of HomingParam(endSwitch, homeSwitch, homeSwitchEdge, indexPulse, direction, hardStop)

endSwitch: float

Do we have an end switch? If so at which end?

homeSwitch: float

Do we have a home switch? If so at which end?

homeSwitchEdge: float

Home switch edge.

indexPulse: bool

Do we have index pulses?

direction: float

Which direction to home to.

hardStop: bool

Perform hard stop homing. End / home switch and index pulse do not have an effect then.

HOMING_METHODS: Dict[being.can.cia_402.HomingParam, int]

CiA 402 homing method lookup.

determine_homing_method(endSwitch: float = 0.0, homeSwitch: float = 0.0, homeSwitchEdge: float = 0.0, indexPulse: bool = False, direction: float = 0.0, hardStop: bool = False) int[source]

Determine homing method number.

Parameters
  • endSwitch (optional) – Do we have an end switch? If so at which end? Default is UNAVAILABLE.

  • homeSwitch (optional) – Do we have a home switch? If so at which end? Default is UNAVAILABLE.

  • homeSwitchEdge (optional) – Home switch edge. Default is UNDEFINED.

  • indexPulse (optional) – Do we have index pulses? Default is False.

  • direction (optional) – Which direction to home to. Default is UNDEFINED.

  • hardStop (optional) – Perform hard stop homing. End / home switch and index pulse do not have an effect then. Default is False.

Returns

Homing method number.

Examples

>>> determine_homing_method()  # Home at current position without moving
35
>>> determine_homing_method(direction=1.0, hardStop=True)  # Forward hard stop homing
-3
>>> determine_homing_method(endSwitch=1.0)  # Forward homing until end switch
18
find_shortest_state_path(start: being.can.cia_402.State, end: being.can.cia_402.State) List[being.can.cia_402.State][source]

Find shortest path from start to end state. Start node is also included in returned path.

Parameters
  • start – Start state.

  • end – Target end state.

Returns

Path from start to end. Empty list for impossible transitions.

Examples

>>> find_shortest_state_path(State.SWITCH_ON_DISABLED, State.OPERATION_ENABLED)
[<State.SWITCH_ON_DISABLED: 3>,
 <State.READY_TO_SWITCH_ON: 4>,
 <State.SWITCHED_ON: 5>,
 <State.OPERATION_ENABLED: 6>]
>>> find_shortest_state_path(State.OPERATION_ENABLED, State.SWITCH_ON_DISABLED)
[<State.OPERATION_ENABLED: 6>, <State.SWITCH_ON_DISABLED: 3>]
>>> find_shortest_state_path(State.OPERATION_ENABLED, State.NOT_READY_TO_SWITCH_ON)
[]  # Not possible to get to NOT_READY_TO_SWITCH_ON!
target_reached(statusword: int) bool[source]

Check if target has been reached from statusword.

Parameters

statusword – Statusword value.

Returns

If target has been reached.

maybe_int(string: str) Union[int, str][source]

Try to cast string to int.

Parameters

string – Input string.

Returns

Maybe an int. Pass on input string otherwise.

Example

>>> maybe_int('123')
123
>>> maybe_int('  0x7b')
123
WHERE_TO_GO_NEXT: Dict[Tuple[being.can.cia_402.State, being.can.cia_402.State], being.can.cia_402.State] = {(<State.START: 1>, <State.NOT_READY_TO_SWITCH_ON: 2>): <State.NOT_READY_TO_SWITCH_ON: 2>, (<State.START: 1>, <State.SWITCH_ON_DISABLED: 3>): <State.NOT_READY_TO_SWITCH_ON: 2>, (<State.START: 1>, <State.READY_TO_SWITCH_ON: 4>): <State.NOT_READY_TO_SWITCH_ON: 2>, (<State.START: 1>, <State.SWITCHED_ON: 5>): <State.NOT_READY_TO_SWITCH_ON: 2>, (<State.START: 1>, <State.OPERATION_ENABLED: 6>): <State.NOT_READY_TO_SWITCH_ON: 2>, (<State.START: 1>, <State.QUICK_STOP_ACTIVE: 7>): <State.NOT_READY_TO_SWITCH_ON: 2>, (<State.NOT_READY_TO_SWITCH_ON: 2>, <State.SWITCH_ON_DISABLED: 3>): <State.SWITCH_ON_DISABLED: 3>, (<State.NOT_READY_TO_SWITCH_ON: 2>, <State.READY_TO_SWITCH_ON: 4>): <State.SWITCH_ON_DISABLED: 3>, (<State.NOT_READY_TO_SWITCH_ON: 2>, <State.SWITCHED_ON: 5>): <State.SWITCH_ON_DISABLED: 3>, (<State.NOT_READY_TO_SWITCH_ON: 2>, <State.OPERATION_ENABLED: 6>): <State.SWITCH_ON_DISABLED: 3>, (<State.NOT_READY_TO_SWITCH_ON: 2>, <State.QUICK_STOP_ACTIVE: 7>): <State.SWITCH_ON_DISABLED: 3>, (<State.SWITCH_ON_DISABLED: 3>, <State.READY_TO_SWITCH_ON: 4>): <State.READY_TO_SWITCH_ON: 4>, (<State.SWITCH_ON_DISABLED: 3>, <State.SWITCHED_ON: 5>): <State.READY_TO_SWITCH_ON: 4>, (<State.SWITCH_ON_DISABLED: 3>, <State.OPERATION_ENABLED: 6>): <State.READY_TO_SWITCH_ON: 4>, (<State.SWITCH_ON_DISABLED: 3>, <State.QUICK_STOP_ACTIVE: 7>): <State.READY_TO_SWITCH_ON: 4>, (<State.READY_TO_SWITCH_ON: 4>, <State.SWITCH_ON_DISABLED: 3>): <State.SWITCH_ON_DISABLED: 3>, (<State.READY_TO_SWITCH_ON: 4>, <State.SWITCHED_ON: 5>): <State.SWITCHED_ON: 5>, (<State.READY_TO_SWITCH_ON: 4>, <State.OPERATION_ENABLED: 6>): <State.SWITCHED_ON: 5>, (<State.READY_TO_SWITCH_ON: 4>, <State.QUICK_STOP_ACTIVE: 7>): <State.SWITCHED_ON: 5>, (<State.SWITCHED_ON: 5>, <State.SWITCH_ON_DISABLED: 3>): <State.SWITCH_ON_DISABLED: 3>, (<State.SWITCHED_ON: 5>, <State.READY_TO_SWITCH_ON: 4>): <State.READY_TO_SWITCH_ON: 4>, (<State.SWITCHED_ON: 5>, <State.OPERATION_ENABLED: 6>): <State.OPERATION_ENABLED: 6>, (<State.SWITCHED_ON: 5>, <State.QUICK_STOP_ACTIVE: 7>): <State.OPERATION_ENABLED: 6>, (<State.OPERATION_ENABLED: 6>, <State.SWITCH_ON_DISABLED: 3>): <State.SWITCH_ON_DISABLED: 3>, (<State.OPERATION_ENABLED: 6>, <State.READY_TO_SWITCH_ON: 4>): <State.READY_TO_SWITCH_ON: 4>, (<State.OPERATION_ENABLED: 6>, <State.SWITCHED_ON: 5>): <State.SWITCHED_ON: 5>, (<State.OPERATION_ENABLED: 6>, <State.QUICK_STOP_ACTIVE: 7>): <State.QUICK_STOP_ACTIVE: 7>, (<State.QUICK_STOP_ACTIVE: 7>, <State.SWITCH_ON_DISABLED: 3>): <State.SWITCH_ON_DISABLED: 3>, (<State.QUICK_STOP_ACTIVE: 7>, <State.READY_TO_SWITCH_ON: 4>): <State.SWITCH_ON_DISABLED: 3>, (<State.QUICK_STOP_ACTIVE: 7>, <State.SWITCHED_ON: 5>): <State.OPERATION_ENABLED: 6>, (<State.QUICK_STOP_ACTIVE: 7>, <State.OPERATION_ENABLED: 6>): <State.OPERATION_ENABLED: 6>, (<State.FAULT_REACTION_ACTIVE: 8>, <State.SWITCH_ON_DISABLED: 3>): <State.FAULT: 9>, (<State.FAULT_REACTION_ACTIVE: 8>, <State.READY_TO_SWITCH_ON: 4>): <State.FAULT: 9>, (<State.FAULT_REACTION_ACTIVE: 8>, <State.SWITCHED_ON: 5>): <State.FAULT: 9>, (<State.FAULT_REACTION_ACTIVE: 8>, <State.OPERATION_ENABLED: 6>): <State.FAULT: 9>, (<State.FAULT_REACTION_ACTIVE: 8>, <State.QUICK_STOP_ACTIVE: 7>): <State.FAULT: 9>, (<State.FAULT_REACTION_ACTIVE: 8>, <State.FAULT: 9>): <State.FAULT: 9>, (<State.FAULT: 9>, <State.SWITCH_ON_DISABLED: 3>): <State.SWITCH_ON_DISABLED: 3>, (<State.FAULT: 9>, <State.READY_TO_SWITCH_ON: 4>): <State.SWITCH_ON_DISABLED: 3>, (<State.FAULT: 9>, <State.SWITCHED_ON: 5>): <State.SWITCH_ON_DISABLED: 3>, (<State.FAULT: 9>, <State.OPERATION_ENABLED: 6>): <State.SWITCH_ON_DISABLED: 3>, (<State.FAULT: 9>, <State.QUICK_STOP_ACTIVE: 7>): <State.SWITCH_ON_DISABLED: 3>}

Lookup for the next intermediate state for a given state transition.

class CiA402Node(nodeId: int, objectDictionary: canopen.objectdictionary.ObjectDictionary, network: canopen.network.Network)[source]

Bases: canopen.node.remote.RemoteNode

Remote CiA 402 node. Communicates with and controls remote drive. Default PDO configuration. State switching helpers. Controlword & statusword communication can happen via SDO or PDO (how argument, 'sdo' and 'pdo').

Caution

Using SDO and PDO for state switching at the same time can lead to problems. E.g. only sending a command via SDO but not setting the same command in the PDO. The outdated PDO value will then interfere when send the next time.

Hint

If the node is constantly in State.NOT_READY_TO_SWITCH_ON, this could indicate deactivated PDO communication. (Default statusword value in PDO is zero which maps to State.NOT_READY_TO_SWITCH_ON).

Note

canopen also has a CiA 402 node implementation (canopen.profiles.p402.BaseNode402). Implemented our own because we wanted more control over SDO / PDO communication and at the time of writing OperationMode.CYCLIC_SYNCHRONOUS_POSITION was not fully supported.

Parameters
  • nodeId – CAN node id to connect to.

  • objectDictionary – Object dictionary for the remote drive.

  • network – Connected network. Mandatory for configuring PDOs during initialization.

setup_txpdo(nr: int, *variables: Union[int, str], overwrite: bool = True, enabled: bool = True, trans_type: being.can.definitions.TransmissionType = TransmissionType.SYNCHRONOUS_CYCLIC, event_timer: Optional[int] = None)[source]

Setup single transmission PDO of node (receiving PDO messages from remote node). Note: Sending / receiving direction always from the remote nodes perspective. Setting event_timer to 0 can lead to KeyErrors on some controllers.

Parameters
  • nr – TxPDO number (1-4).

  • *variables – CANopen variables to register to receive from remote node via TxPDO.

  • enabled – Enable or disable TxPDO.

  • overwrite – Overwrite TxPDO.

  • trans_type – Event based or synchronized transmission

  • event_timer

setup_rxpdo(nr: int, *variables: Union[int, str], overwrite: bool = True, enabled: bool = True, trans_type: being.can.definitions.TransmissionType = TransmissionType.SYNCHRONOUS_CYCLIC)[source]

Setup single receiving PDO of node (sending PDO messages to remote node). Note: Sending / receiving direction always from the remote nodes perspective.

Parameters
  • nr – RxPDO number (1-4).

  • *variables – CANopen variables to register to send to remote node via RxPDO.

  • enabled – Enable or disable RxPDO.

  • overwrite – Overwrite RxPDO.

  • trans_type – Event based or synchronized transmission

get_state(how: str = 'sdo') being.can.cia_402.State[source]

Get current node state.

Parameters

how (optional) – Which communication channel to use. Either via 'sdo' or 'pdo'. 'sdo' by default.

Returns

Current CiA 402 state.

set_state(target: being.can.cia_402.State, how: str = 'sdo')[source]

Set node to a new target state. Target state has to be reachable from node’s current state. RuntimeError otherwise.

Parameters
  • target – Target state to switch to.

  • how (optional) – Communication channel. 'sdo' (default) or 'pdo'.

state_switching_job(target: being.can.cia_402.State, how: str = 'sdo', timeout: float = 1.0) Iterator[being.can.cia_402.State][source]

Create a state switching job generator. The generator will check the current state during each cycle and steer the state machine towards the desired target state (traversing necessary intermediate accordingly). Implemented as generator so that multiple nodes can be switched in parallel.

Parameters
  • target – Target state to switch to.

  • how (optional) – Communication channel. 'sdo' (default) or 'pdo'.

  • timeout (optional) – Optional timeout value in seconds. 1.0 second by default.

Yields

Current states.

change_state(target: being.can.cia_402.State, how: str = 'sdo', timeout: float = 1.0) Union[being.can.cia_402.State, Iterator[being.can.cia_402.State]][source]

Change to a specific target state and traverse necessary intermediate states. Blocking.

Parameters
  • target – Target state to switch to.

  • how (optional) – Communication channel. 'sdo' (default) or 'pdo'.

  • timeout (optional) – Optional timeout value in seconds. 1.0 second by default.

Returns

Final state.

get_operation_mode() being.can.cia_402.OperationMode[source]

Get current operation mode.

set_operation_mode(op: being.can.cia_402.OperationMode)[source]

Set operation mode.

Parameters

op – New target mode of operation.

restore_states_and_operation_mode(how='sdo', timeout: float = 2.0)[source]

Restore NMT state, CiA 402 state and operation mode. Implemented as context manager.

Parameters
  • how (optional) – Communication channel. 'sdo' (default) or 'pdo'.

  • timeout (optional) – Timeout duration.

Example

>>> with node.restore_states_and_operation_mode():
...     # Do something fancy with the states
...     pass

Warning

Deprecated. Led to more problems than it solved…

reset_fault()[source]

Perform fault reset to SWITCH_ON_DISABLED.

switch_off(timeout: float = 1.0)[source]

Switch off drive. Same state as on power-up.

Parameters

timeout (optional) – Timeout duration.

disable(timeout: float = 1.0)[source]

Disable drive (no power).

Parameters

timeout (optional) – Timeout duration.

enable(timeout: float = 1.0)[source]

Enable drive.

Parameters

timeout (optional) – Timeout duration.

set_target_position(pos)[source]

Set target position in device units.

get_actual_position()[source]

Get actual position in device units.

set_target_velocity(vel)[source]

Set target velocity in device units.

get_actual_velocity()[source]

Get actual velocity in device units.

move_to(position: int, velocity: Optional[int] = None, acceleration: Optional[int] = None, immediately: bool = True)[source]

Move to position. For OperationMode.PROFILED_POSITION.

Parameters
  • position – Target position.

  • velocity – Profile velocity (if any).

  • acceleration – Profile acceleration / deceleration (if any).

  • immediately – If True overwrite ongoing command.

move_with(velocity: int, acceleration: Optional[int] = None, immediately: bool = True)[source]

Move with velocity. For OperationMode.PROFILE_VELOCITY.

Parameters
  • velocity – Target velocity.

  • acceleration – Profile acceleration / deceleration (if any).

  • immediately – If True overwrite ongoing command.

manufacturer_device_name()[source]

Get manufacturer device name.

apply_settings(settings: Dict[str, Any])[source]

Apply multiple settings to CANopen node. Path syntax for nested entries but it is also possible to use numbers, bin and hex notation for path entries. E.g. someName/0x00 (see maybe_int()).

Parameters

settings – Settings to apply. Addresses (path syntax) -> value entries.

Example

>>> settings = {
...     'Software Position Limit/Minimum Position Limit': 0,
...     'Software Position Limit/Maximum Position Limit': 10000,
... }
... node.apply_settings(settings)

being.can.definitions module

Some CANopen definitions.

class FunctionCode(value)[source]

Bases: enum.IntEnum

Canopen function operation codes.

Todo

Is FunctionCode the right name for this?

NMT = 0x0

0x0 + node id

SYNC = 0x80

0x80 + node id

EMERGENCY = 0x80

0x80 + node id

PDO1tx = 0x180

0x180 + node id

PDO1rx = 0x200

0x200 + node id

PDO2tx = 0x280

0x280 + node id

PDO2rx = 0x300

0x300 + node id

PDO3tx = 0x380

0x380 + node id

PDO3rx = 0x400

0x400 + node id

PDO4tx = 0x480

0x480 + node id

PDO4rx = 0x500

0x500 + node id

SDOtx = 0x580

0x580 + node id

SDOrx = 0x600

0x600 + node id

NMTErrorControl = 0x700

0x700 + node id

class TransmissionType(value)[source]

Bases: enum.IntEnum

PDO transmission type.

SYNCHRONOUS_ACYCLIC = 0
SYNCHRONOUS_CYCLIC = 1
SYNCHRONOUS_RTR = 252
ASYNCHRONOUS_RTR = 253
ASYNCHRONOUS_INTERNAL = 254
ASYNCHRONOUS = 255

being.can.nmt module

NMT states. String constants for the canopen NMT commands.

OPERATIONAL: str = 'OPERATIONAL'

All CANopen services can be used.

STOPPED: str = 'STOPPED'

No CANopen services can be used, except NMT and Heartbeat.

SLEEP: str = 'SLEEP'

Newer CiA 320 NMT state?

PRE_OPERATIONAL: str = 'PRE-OPERATIONAL'

All CANopen services can be used, except PDO services.

INITIALISING: str = 'INITIALISING'

Node is initialising.

RESET: str = 'RESET'

Reset.

RESET_COMMUNICATION: str = 'RESET COMMUNICATION'

Reset communication. Can be used to resolve PDO communication errors.

being.can.pcan_darwin_patch module

Temporary workaround for a small bug when using python-can on a Mac with a PCAN interface running with libPCBUSB == 0.9. More details can be found here: https://github.com/hardbyte/python-can/issues/957.

Caution

This issue seems to be fixed with python-can version >= 4.0.0. See https://github.com/hardbyte/python-can/blob/develop/CHANGELOG.md

is_pcan_lib_installed() bool[source]

Check if PCAN driver library is installed or not.

does_python_can_need_patching() bool[source]

Check python-can version number for issue.

patch_pcan_on_darwin()[source]

Temporary workaround for an issue with the PCAN interface on a Mac and libPCBUSB version 0.9 (32/64 bit data type issue). Patches PCAN message structures in python-can (can.interfaces.pcan).

Example

>>> import can
... import canopen
... # Import can & canopen before patching
... patch_pcan_on_darwin()